Skip to content

Conversation

@Pitrified
Copy link

Thanks to https://answers.gazebosim.org/question/12118/intermittent-segmentation-fault-possibly-by-custom-worldplugin-attaching-and-detaching-child/?answer=24271#post-id-24271

If the call to Detach is done during an update of the physics engine, a
joint that was present in the beginning of the iteration of the physics
engine is suddenly erased by the call to the Detach function, resulting
in a segmentation fault.

The solution is to save the joints in a vector during the detach_callback,
and execute the actual Detach in another callback, linked to the event
ConnectBeforePhysicsUpdate.

Thanks to https://answers.gazebosim.org/question/12118/intermittent-segmentation-fault-possibly-by-custom-worldplugin-attaching-and-detaching-child/?answer=24271#post-id-24271

If the call to Detach is done during an update of the physics engine, a
joint that was present in the beginning of the iteration of the physics
engine is suddenly erased by the call to the Detach function, resulting
in a segmentation fault.

The solution is to save the joints in a vector during the detach_callback,
and execute the actual Detach in another callback, linked to the event
ConnectBeforePhysicsUpdate.
@awesomebytes
Copy link
Collaborator

awesomebytes commented Apr 29, 2020

That's a great contribution, thanks @Pitrified!

I did experience some isolated random crashes some times and I had no clue why, this makes a lot of sense.

I don't have time to try it right now, but I'll give it a try and merge it when I do (in a month maybe).

@idoria75
Copy link

idoria75 commented May 3, 2020

I can recommend the solution provided by @Pitrified. I have been using the plugin almost every day for the last 6 months and my simulation would crash quite often as I perform multiple detaches in different times during my scenario. The crashes were gone after applying the solution provided by bwibrin (4 months of daily usage now).

One thing to note: The crashes may happen again if Island Threads are being used, though not as often as before. Haven't found a solution for this yet, but will update here if I find a solution for that.

@awesomebytes
Copy link
Collaborator

@idoria75 thanks for the great feedback. I still need a bit of time to build, run and play around with it at some point. I actually would like to be to reproduce the bug automatically somehow (stressing a lot a simple example?) and then see how it doesn't happen anymore after this patch (which I totally believe it works).

@idoria75
Copy link

idoria75 commented May 3, 2020

@awesomebytes of course, take your time. I just wanted to share my experience using the plugin and also mention the issue with multithreading. I spent a couple of weeks trying to figure out the issue/fix myself but could never really fix it before the mentioned solution came up.

Unfortunately I don't have my test case to share anymore, but if you would like a hand on that, I could try to replicate a similar situation using the provided demo scenario. As it has been of great use to me, it's only fair that I can offer something back somehow.

@Dale-Koenig
Copy link

Worked for me. Spamming detach/attach, it would crash maybe one in 20-30 times before, and hasn't crashed since this fix.

Comment on lines +18 to +19
std::vector<fixedJoint> vect;
this->detach_vector = vect;
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't think this is necessary.

fixedJoint j;
if(this->getJoint(model1, link1, model2, link2, j)){
j.joint->Detach();
this->detach_vector.push_back(j);
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I believe this operation should be protected by a mutex.

If I understand correctly, the cause of the crash is that sometimes the detach operation was called during the physics update loop, that's why you must postpone it and do it in later in the update callback.

Then it is possible that you are both reading and writing on the vector at the same time, and should be protected by a mutex.

// thanks to https://answers.gazebosim.org/question/12118/intermittent-segmentation-fault-possibly-by-custom-worldplugin-attaching-and-detaching-child/?answer=24271#post-id-24271
void GazeboRosLinkAttacher::OnUpdate()
{
if(!this->detach_vector.empty())
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This should also be protected by a mutex for the reason above.

guptavaibhav0 added a commit to epfl-lasa/gazebo_ros_link_attacher that referenced this pull request Dec 17, 2020
yizhengzhang1 pushed a commit to yizhengzhang1/gazebo_ros_link_attacher that referenced this pull request Aug 21, 2021
yizhengzhang1 pushed a commit to yizhengzhang1/gazebo_ros_link_attacher that referenced this pull request Aug 21, 2021
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

5 participants